Skip to content

QOS Profile support#1150

Open
Roald-Schaum wants to merge 13 commits intoRobotWebTools:ros2from
SHC-ASTRA:ros2
Open

QOS Profile support#1150
Roald-Schaum wants to merge 13 commits intoRobotWebTools:ros2from
SHC-ASTRA:ros2

Conversation

@Roald-Schaum
Copy link

@Roald-Schaum Roald-Schaum commented Feb 18, 2026

Public API Changes

register_advertisement now has a QoSProfile variable named 'qos'
subscribe now has a QoSProfile variable named 'qos'

If the qos variable is not supplied at any point in the pipeline, it defaults to the currently preexisting QOS settings.

Description

Message topics now have support for QOS profiles. This was not a thing in ROS1, but with ROS 2 it is necessary to have compliant QOS profiles between all publishers and subscribers on a node.

#887

@Roald-Schaum Roald-Schaum marked this pull request as draft February 18, 2026 02:35
@Roald-Schaum Roald-Schaum marked this pull request as ready for review February 18, 2026 03:50
@bjsowa
Copy link
Member

bjsowa commented Mar 4, 2026

Thank you for the PR! QoS support has been a long awaited feature in Rosbridge. As this is extending the protocol, it will need more thorough discussion on the changes. I summon @EzraBrooks @MatthijsBurgh @sea-bass .

In the meantime, could you update the Protocol Specification file (ROSBRIDGE_PROTOCOL.md) ?

@Roald-Schaum
Copy link
Author

I sincerely apologize for how many commits this has been, I can't actually test any of the code on my own system because of a very abnormal ROS setup that I have, so I've been relying on the github actions to verify if my code actually works.

@Roald-Schaum
Copy link
Author

These tests failures are from the tests having incompatible QoS settings between the publishers and subscribers. They all pass if the change is made, but wasn't sure if it is my place to change them.

@MatthijsBurgh
Copy link
Contributor

I have seen this PR. I will try to review as soon as possible. But probably require 1 week.

Comment on lines +223 to +231
# Shouldn't need to attempt this now
# infos = self.node_handle.get_publishers_info_by_topic(self.topic)

# if len(infos) > 0 and all(
# pub.qos_profile.durability == DurabilityPolicy.TRANSIENT_LOCAL for pub in infos
# ):
# self.qos.durability = DurabilityPolicy.TRANSIENT_LOCAL
# if any(pub.qos_profile.reliability == ReliabilityPolicy.BEST_EFFORT for pub in infos):
# self.qos.reliability = ReliabilityPolicy.BEST_EFFORT
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

remove commented code

Comment on lines +381 to +382
* **qos** - the qos profile of the topic to subscribe to. If not specified,
queue_depth is set to 10
Copy link
Contributor

@EzraBrooks EzraBrooks Mar 5, 2026

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

If we're already changing the default queue depth from 100 to 10, I would argue we should break the convention entirely and use a QoSProfile object (defaulting to the default QoS) for this state internally instead of that strange QoSProfile | int type.

Copy link
Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I agree that it's strange, but that's what the official rclpy docs use.

The reason I changed the default queue_depth to 10 is because of the QoS wiki entry kilted (also on rolling) states that is the default queue_depth. I'm open to changing those back, and removing the QoSProfile | int type, but I figured I'd try to make it more consistent with the more easily accessed docs.

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I'm more concerned about the strange union type than I am about the change in the default value, to be honest

(optional) "fragment_size": <int>,
(optional) "compression": <string>
(optional) "compression": <string>,
(optional) "qos": <QoSProfile>
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This doesn't really correspond to how the qos is retrieved in the implementation, where you try to resolve the qos_depth, durability_policy, etc.

Though, IMO it would look better as a nested structure, for example qos.depth, qos.durability, etc.

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment

Labels

None yet

Projects

None yet

Development

Successfully merging this pull request may close these issues.

4 participants